roscpp overview: Initialization and Shutdown | Basics | Advanced: Traits [ROS C Turtle] | Advanced: Custom Allocators [ROS C Turtle] | Advanced: Serialization and Adapting Types [ROS C Turtle] | Publishers and Subscribers | Services | Parameter Server | Timers (Periodic Callbacks) | NodeHandles | Callbacks and Spinning | Logging | Names and Node Information | Time | Exceptions | Compilation Options | Advanced: Internals | tf/Overview | tf/Tutorials | C++ Style Guide

roscpp 不会去尝试为你的应用指定一个线程模型。这意味着尽管roscpp可能会在后台使用线程进行网络管理、安排调度或者其他一些工作,它也始终不会将自己的线程暴露给你的应用(就是说它是不会让你用它的线程进行用户定义的工作的)。但是,如果你愿意,roscpp允许你的回调函数从任意数量的线程中被调用。接下来的教程将会指导你开设线程,并在线程中开始调用你的回调函数。

最终的结果是你需要进行一些线程调度与配置工作,才能让你的订阅、你的服务或者其他的回调工作能够被正确的调用。最常用的解决方案是使用 ros::spin(), 不过你也可以选择使用下述的其他选项之一。

注意: 回调的队列/轮询不会对roscpp内部的网络通信产生任何影响。它们只会在用户的回调发生时产生作用。它们将会对订阅队列产生一个影响,这个影响取决于你处理回调的速度以及消息到来的速度,这些速度的快慢将会决定是否有消息会被丢弃。

单线程轮询

首先我们考虑一种最简单也最为常用的情况,最简单也最为常用的单线程轮询方式是使用ros::spin()

   1 ros::init(argc, argv, "my_node");
   2 ros::NodeHandle nh;
   3 ros::Subscriber sub = nh.subscribe(...);
   4 ...
   5 ros::spin();

在这个简单的应用中,所有的用户回调都会在ros::spin()内部被调用。 ros::spin() 将会一直工作直到它所在的节点被关闭,关闭的方式有调用ros::shutdown() 或者在终端按下 Ctrl-C.

另一种常见的方式是周期性地调用 ros::spinOnce()

   1 ros::Rate r(10); // 10 hz
   2 while (should_continue)
   3 {
   4   ... do some work, publish some messages, etc. ...
   5   ros::spinOnce();
   6   r.sleep();
   7 }

ros::spinOnce() 将会在某一个时间点上调用所有正在等待中的回调函数。

当然,我们自己也是可以来实现一个spin()的,这个也很简单,参考下面的代码:

   1 #include <ros/callback_queue.h>
   2 ros::NodeHandle n;
   3 while (ros::ok())
   4 {
   5   ros::getGlobalCallbackQueue()->callAvailable(ros::WallDuration(0.1));
   6 }

上面这个代码的意思是:以0.1秒的时间间隔进行轮询,等待回调函数被调用。

编写一个自己的spinOnce()也很简单,只要将ros::WallDuration()中的时间间隔设置为0即可:

   1 #include <ros/callback_queue.h>
   2 
   3 ros::getGlobalCallbackQueue()->callAvailable(ros::WallDuration(0));

注意: spin()spinOnce()是为单线程应用而设计的,在多线程的调用中没有被优化。如果你的应用中需要在多线程中进行轮询,那么请看下面的多线程轮询章节。

多线程轮询

roscpp provides some built-in support for calling callbacks from multiple threads. There are two built-in options for this:

ros::MultiThreadedSpinner

  • MultiThreadedSpinner is a blocking spinner, similar to ros::spin(). You can specify a number of threads in its constructor, but if unspecified (or set to 0), it will use a thread for each CPU core.

       1 ros::MultiThreadedSpinner spinner(4); // Use 4 threads
       2 spinner.spin(); // spin() will not return until the node has been shutdown
       3 
    

ros::AsyncSpinner (since 0.10)

  • AsyncSpinner API (Jade)

  • A more useful threaded spinner is the AsyncSpinner. Instead of a blocking spin() call, it has start() and stop() calls, and will automatically stop when it is destroyed. An equivalent use of AsyncSpinner to the MultiThreadedSpinner example above, is:

       1 ros::AsyncSpinner spinner(4); // Use 4 threads
       2 spinner.start();
       3 ros::waitForShutdown();
    
  • Please note that the ros::waitForShutdown() function does not spin on its own, so the example above will spin with 4 threads in total.

CallbackQueue::callAvailable() and callOne()

See also: CallbackQueue API docs

You can create callback queues this way:

#include <ros/callback_queue.h>
...
ros::CallbackQueue my_queue;

The CallbackQueue class has two ways of invoking the callbacks inside it: callAvailable() and callOne(). callAvailable() will take everything currently in the queue and invoke all of them. callOne() will simply invoke the oldest callback on the queue.

Both callAvailable() and callOne() can take in an optional timeout, which is the amount of time they will wait for a callback to become available before returning. If this is zero and there are no callbacks in the queue the method will return immediately.

Through ROS 0.10 the default timeout has been 0.1 seconds. ROS 0.11 makes the default 0.

Advanced: Using Different Callback Queues

You may have noticed the call to ros::getGlobalCallbackQueue() in the above implementation of spin(). By default, all callbacks get assigned into that global queue, which is then processed by ros::spin() or one of the alternatives. roscpp also lets you assign custom callback queues and service them separately. This can be done in one of two granularities:

  1. Per subscribe(), advertise(), advertiseService(), etc.

  2. Per NodeHandle

(1) is possible using the advanced versions of those calls that take a *Options structure. See the API docs for those calls for more information.

(2) is the more common way:

   1 ros::NodeHandle nh;
   2 nh.setCallbackQueue(&my_callback_queue);

This makes all subscription, service, timer, etc. callbacks go through my_callback_queue instead of roscpp's default queue. This means ros::spin() and ros::spinOnce() will not call these callbacks. Instead, you must service that queue separately. You can do so manually using the ros::CallbackQueue::callAvailable() and ros::CallbackQueue::callOne() methods:

   1 my_callback_queue.callAvailable(ros::WallDuration());
   2 // alternatively, .callOne(ros::WallDuration()) to only call a single callback instead of all available
   3 

The various *Spinner objects can also take a pointer to a callback queue to use rather than the default one:

   1 ros::AsyncSpinner spinner(0, &my_callback_queue);
   2 spinner.start();

or

   1 ros::MultiThreadedSpinner spinner(0);
   2 spinner.spin(&my_callback_queue);

Uses

Separating out callbacks into different queues can be useful for a number of reasons. Some examples include:

  1. Long-running services. Assigning a service its own callback queue that gets serviced in a separate thread means that service is guaranteed not to block other callbacks.
  2. Threading specific computationally expensive callbacks. Similar to the long-running service case, this allows you to thread specific callbacks while keeping the simplicity of single-threaded callbacks for the rest your application.

    ——翻译工作尚未结束,我会在后续陆续完成本章的翻译工作。也希望更多的ros爱好者加入翻译工作中,用我们的双手去创造中国机器人事业的未来:github id: HaskiDuan——

Wiki: roscpp/Overview/Callbacks and Spinning/cn (last edited 2017-08-26 11:48:32 by huskyduan)